Digital Twin Troubleshooting
Physics parameters
Object slipping from multi-finger gripper
Problem: I have a robot configured with a mutli-finger gripper, but after closing the gripper and moving the arm, the object slips from its fingers.
Solution: Increase impratio
and enable multiccd
for more information read Preventing slip:
<option integrator="implicitfast">
<flag multiccd="enable" />
</option>
<option cone="elliptic" impratio="10" />
Error: mass and inertia of moving bodies must be larger than mjMINVAL
Problem: When launching MoveIt Pro, it fails to launch with an error message "mass and inertia of moving bodies must be larger than mjMINVAL".
The following example is a link missing inertial values
WARNING: Geom with duplicate name '' encountered in URDF, creating an unnamed geom.
Error: mass and inertia of moving bodies must be larger than mjMINVAL
Element name 'wrist_link', id 11
The warning can be ignored, and the issue with mjMINVAL is because the link does not specify any inertia, which mujoco interprets as 0.
Solution: Add inertial values:
Change
<link name="wrist_link"/>
To
<link name="wrist_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.05"/>
<inertia ixx="1.0E-05" ixy="0" ixz="0" iyy="1.0E-05" iyz="0" izz="1.0E-05"/>
</inertial>
</link>
Robot arm struggles to achieve expected movement
Problem: When I command motion for my robot, the movement is slow or weak and may not achieve the goal.
Solution: If the robot is very weak, incorrect actuator force limits may have been set in the urdf.
This can happen if the URDF uses different units or scale than MJCF.
Remove “actuatorfrcrange” statements from XML - these limit the actuator force range actuatorfrcrange="-20 20"
.
Robot arm is jittery and unable to move
Problem: When the robot is idle or being commanded a motion, the robot is jittery and unable to move.
Solution: Your actuator Kp may be too high, and the simulation is resetting. Try adjusting the following values:
<position
class="robot"
name="linear_rail_joint"
joint="linear_rail_joint"
kp="750"
dampratio="1.0"
/>
Robot description
Xacro arguments are not parsed properly
Problem: Xacro arguments are not parsed properly.
Solution: Refer to our Xacro Troubleshooting page here.
Error: number of faces should be between 1 and 200000
Problem: When launching MoveIt Pro, it fails to launch with an error message involving "number of faces".
Error: number of faces should be between 1 and 200000 in STL file '../../body.stl'; perhaps this is an ASCII file?
Element name 'body', id 0
Solution: You may need to git lfs pull
, but if the STL file actually does have more than 200,000 faces, you can reduce the number of faces (the resolution of the object) in the STL file using the following script decimate.sh
:
./decimate.sh body.stl body_decimated.stl
#!/bin/bash
# decimate_mesh.sh
# A Bash script to decimate an STL mesh to 10% of its original face count using Blender.
# Exit immediately if a command exits with a non-zero status.
set -e
# Function to display usage information
usage() {
echo "Usage: $0 input_file.stl output_file.stl"
echo "Example: $0 model_original.stl model_decimated.stl"
exit 1
}
# Check if exactly two arguments are provided
if [ "$#" -ne 2 ]; then
echo "Error: Incorrect number of arguments."
usage
fi
# Assign input and output file paths
INPUT_FILE="$1"
OUTPUT_FILE="$2"
# Check if input file exists
if [ ! -f "$INPUT_FILE" ]; then
echo "Error: Input file '$INPUT_FILE' does not exist."
exit 1
fi
# Check if Blender is installed
if ! command -v blender &> /dev/null; then
echo "Error: Blender is not installed or not found in PATH."
exit 1
fi
# Inform the user that the decimation process is starting
echo "Decimating '$INPUT_FILE' to '$OUTPUT_FILE' with 10% of the original faces..."
# Execute Blender in background mode with an embedded Python script
blender --background --python-exit-code 1 --python /dev/stdin -- "$INPUT_FILE" "$OUTPUT_FILE" <<EOF
import bpy
import sys
def main():
# Retrieve input and output file paths from command-line arguments
argv = sys.argv
if "--" not in argv:
print("Usage: blender --background --python script.py -- input.stl output.stl")
sys.exit(1)
idx = argv.index("--")
if len(argv) < idx + 3:
print("Error: Not enough arguments provided.")
sys.exit(1)
input_file = argv[idx + 1]
output_file = argv[idx + 2]
# Clear existing objects
bpy.ops.wm.read_factory_settings(use_empty=True)
# Import the STL file
bpy.ops.import_mesh.stl(filepath=input_file)
# Assume the imported object is the active object
obj = bpy.context.selected_objects[0]
bpy.context.view_layer.objects.active = obj
# Switch to Object Mode
bpy.ops.object.mode_set(mode='OBJECT')
# Apply the Decimate modifier
decimate_modifier = obj.modifiers.new(name="Decimate", type='DECIMATE')
decimate_modifier.ratio = 0.10 # Reduce to 10% of original faces
decimate_modifier.use_collapse_triangulate = True # Optional: Triangulate after decimation
# Apply the modifier
bpy.ops.object.modifier_apply(modifier=decimate_modifier.name)
# Optional: Recalculate normals to fix any issues
bpy.ops.object.mode_set(mode='EDIT')
bpy.ops.mesh.select_all(action='SELECT')
bpy.ops.mesh.normals_make_consistent(inside=False)
bpy.ops.object.mode_set(mode='OBJECT')
# Export the decimated mesh as STL
bpy.ops.export_mesh.stl(filepath=output_file, use_selection=True)
print(f"Decimation complete. Output saved to '{output_file}'.")
if __name__ == "__main__":
main()
EOF
# Check if Blender executed successfully
if [ "$?" -ne 0 ]; then
echo "Error: Blender encountered an issue during decimation."
exit 1
fi
# Inform the user that the process was successful
echo "Successfully decimated '$INPUT_FILE' to '$OUTPUT_FILE'."
exit 0
After generating the file, find and replace body.stl with body_decimated.stl in all XML files
ros2_control node terminates with "Wrong state or command interface configuration" error
Problem: When launching MoveIt Pro, it fails to launch with an error message involving state or command interfaces.
drivers-1 | [ros2_control_node-1] terminate called after throwing an instance of 'std::runtime_error'
drivers-1 | [ros2_control_node-1] what(): Wrong state or command interface configuration.
drivers-1 | [ros2_control_node-1] missing state interfaces:
drivers-1 | [ros2_control_node-1]
drivers-1 | [ros2_control_node-1] missing command interfaces:
drivers-1 | [ros2_control_node-1] ' yumi_joint_1_l/position ' ' yumi_joint_1_l/velocity ' ' yumi_joint_2_l/position ' ' yumi_joint_2_l/velocity ' ' yumi_joint_7_l/position ' ' yumi_joint_7_l/velocity ' ' yumi_joint_3_l/position ' ' yumi_joint_3_l/velocity '' yumi_joint_4_l/position ' ' yumi_joint_4_l/velocity ' ' yumi_joint_5_l/position ' ' yumi_joint_5_l/velocity ' ' yumi_joint_6_l/position ' ' yumi_joint_6_l/velocity ' ' yumi_joint_1_r/position ' ' yumi_joint_1_r/velocity ' ' yumi_joint_2_r/position ' ' yumi_joint_2_r/velocity ' ' yumi_joint_7_r/position ' ' yumi_joint_7_r/velocity ' ' yumi_joint_3_r/position ' ' yumi_joint_3_r/velocity ' ' yumi_joint_4_r/position ' ' yumi_joint_4_r/velocity ' ' yumi_joint_5_r/position ' ' yumi_joint_5_r/velocity ' ' yumi_joint_6_r/position ' ' yumi_joint_6_r/velocity ' ' gripper_l_joint/position ' ' gripper_l_joint/velocity ' ' gripper_r_joint/position ' ' gripper_r_joint/velocity '
Solution: The mujoco sim sim only simulates velocity or position command interfaces, you cannot create both, which MoveIt Stup Assistant (MSA) does by default. Remove the velocity command_interface from ros_controllers.yaml and your robot's ros2_control xacro:
left_arm_controller:
ros_parameters:
joints:
- yumi_joint_1_l
- yumi_joint_2_l
- yumi_joint_7_l
- yumi_joint_3_l
- yumi_joint_4_l
- yumi_joint_5_l
- yumi_joint_6_l
command_interfaces:
- position
**- velocity**
state_interfaces:
- position
- velocity
allow_nonzero_velocity_at_trajectory_end: true
<joint name="yumi_joint_1_l">
<command_interface name="position"/>
<command_interface name="velocity"/>
<state_interface name="position">
<param name="initial_value">${initial_positions['yumi_joint_1_l']}</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>